Class KeyFrame

Class Documentation

class KeyFrame

Class to store the necessary information of a keyframe, including index, current pose, key points and corresponding descriptors, etc.

Public Functions

KeyFrame() = default
KeyFrame(double _time_stamp, int _index, Vector3d &_vio_T_w_i, Matrix3d &_vio_R_w_i, cv::Mat &_image, vector<cv::Point3f> &_point_3d, vector<cv::Point2f> &_point_2d_uv, vector<cv::Point2f> &_point_2d_normal, vector<double> &_point_id, int _sequence)

New keyframe creation from scratch.

Parameters
  • _time_stamp – New keyframe time stamp.

  • _index – New keyframe index.

  • _vio_T_w_i – New keyframe translation (vector3d) from current pose to global frame.

  • _vio_R_w_i – New keyframe rotation (matrix3d) from current pose to global frame.

  • _image – New keyframe image (for descriptor extraction, released soon).

  • _point_3d – vector of all the 3D key points belonging to this keyframe.

  • _point_2d_uv – vector of all the raw 2D key points belonging to this keyframe.

  • _point_2d_normal – vector of all the homogeneous undistorted 2D key points belonging to this keyframe.

  • _point_id – vector of the corresponding index of the points.

  • _sequence – current sequence that the new keyframe should belong to.

KeyFrame(double _time_stamp, int _index, Vector3d &_vio_T_w_i, Matrix3d &_vio_R_w_i, Vector3d &_T_w_i, Matrix3d &_R_w_i, cv::Mat &_image, int _loop_index, Eigen::Matrix<double, 8, 1> &_loop_info, vector<cv::KeyPoint> &_keypoints, vector<cv::KeyPoint> &_keypoints_norm, vector<BRIEF::bitset> &_brief_descriptors)

Loaded keyframe from prior pose graph map.

Parameters
  • _time_stamp – Loaded keyframe time stamp.

  • _index – Loaded keyframe index.

  • _vio_T_w_i – Loaded keyframe translation (vector3d) from its pose to initial frame.

  • _vio_R_w_i – Loaded keyframe rotation (matrix3d) from its pose to initial frame.

  • _T_w_i – Loaded keyframe translation (vector3d) from its pose to global frame.

  • _R_w_i – Loaded keyframe rotation (matrix3d) from its pose to global frame.

  • _image – Loaded keyframe image (for descriptor extraction, released soon).

  • _loop_index – The index of its associated old key frame index.

  • _loop_info – The relative transform between current and associated old key frame.

  • _keypoints – Vector of raw key points.

  • _keypoints_norm – Vector of 2D undistorted key points.

  • _brief_descriptors – Vector of corresponding brief descriptors of the key points.

bool findConnection(std::shared_ptr<KeyFrame> &old_kf)

Find the connection thus acquire relative transform between current frame and the loop frame.

Parameters

old_kf – The old keyframe that was detected by PoseGraph::detectLoop.

Returns

True if loop has been detected.

void computeWindowBRIEFPoint()

Compute windowed brief descriptors according to the corresponding key points.

void computeBRIEFPoint()

Compute fast corner detector and corresponding brief descriptors.

int HammingDis(const BRIEF::bitset &a, const BRIEF::bitset &b)

Hamming distance between two BRIEF descriptors to get the similarity.

Returns

Hamming distance.

bool searchInArea(const BRIEF::bitset window_descriptor, const std::vector<BRIEF::bitset> &descriptors_old, const std::vector<cv::KeyPoint> &keypoints_old, const std::vector<cv::KeyPoint> &keypoints_old_norm, cv::Point2f &best_match, cv::Point2f &best_match_norm)

Search the best match index and point given vector of all previous descriptors.

Parameters
  • window_descriptor – Descriptor in a window of the inquiry keyframe.

  • descriptors_old – The vector of old descriptors.

  • keypoints_old – The vector of old keypoints (raw).

  • keypoints_old_norm – The vector of old keypoints (undistorted).

  • best_match[out] Assign the best matched point from keypoints_old.

  • best_match_norm[out] Assign the best matched point from keypoints_old_norm.

Returns

true if a best match has been found; false otherwise.

void searchByBRIEFDes(std::vector<cv::Point2f> &matched_2d_old, std::vector<cv::Point2f> &matched_2d_old_norm, std::vector<uchar> &status, const std::vector<BRIEF::bitset> &descriptors_old, const std::vector<cv::KeyPoint> &keypoints_old, const std::vector<cv::KeyPoint> &keypoints_old_norm)

Generate the collection of best matches according to current and previous 2D points with descriptors.

Parameters
  • matched_2d_old[out] Collection of points belonging to old frames that best match current frame.

  • matched_2d_old_norm[out] Collection of undistorted points belonging to old frames that best match current frame.

  • status[out] Vector of flags representing whether a best match has been found for each point.

  • descriptors_old – The vector of old descriptors, waiting to be compared.

  • keypoints_old – The vector of old keypoints (raw).

  • keypoints_old_norm – The vector of old keypoints (undistorted).

void FundmantalMatrixRANSAC(const std::vector<cv::Point2f> &matched_2d_cur_norm, const std::vector<cv::Point2f> &matched_2d_old_norm, vector<uchar> &status)
void PnPRANSAC(const vector<cv::Point2f> &matched_2d_old_norm, const std::vector<cv::Point3f> &matched_3d, std::vector<uchar> &status, Eigen::Vector3d &PnP_T_old, Eigen::Matrix3d &PnP_R_old)

Get the inliers and pose of old frame features (to be matched).

Parameters
  • matched_2d_old_norm – Vector of 2D image points in image plane.

  • matched_3d – Vector of 3D landmark points in camera coordinate space.

  • status[out] Output vector that represents whether a point is inlier via RANSAC.

  • PnP_T_old[out] Translation vector from old landmark frame to initial frame.

  • PnP_R_old[out] Rotation matrix from old landmark frame to initial frame.

void getVioPose(Eigen::Vector3d &_T_w_i, Eigen::Matrix3d &_R_w_i)

Get the VIO pose of this keyframe.

Parameters
  • _T_w_i[out] Translation vector3d from current vio pose to world.

  • _R_w_i[out] Rotational matrix3d from current vio pose to world.

void getPose(Eigen::Vector3d &_T_w_i, Eigen::Matrix3d &_R_w_i)

Get the pose of this keyframe.

Parameters
  • _T_w_i[out] Translation vector3d from current pose to world.

  • _R_w_i[out] Rotational matrix3d from current pose to world.

void updatePose(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i)

Update pose of the keyframe.

Parameters
  • _T_w_i – Input translation vector3d from current pose to world.

  • _R_w_i – Input rotational matrix3d from current pose to world.

void updatePose_noz(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i)

Update pose of the keyframe ignoring z axis.

Parameters
  • _T_w_i – Input translation vector3d from current pose to world.

  • _R_w_i – Input rotational matrix3d from current pose to world.

void updateVioPose(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i)

Update pose together with VIO pose of the keyframe.

Parameters
  • _T_w_i – Input translation vector3d from current pose to world.

  • _R_w_i – Input rotational matrix3d from current pose to world.

void updateVioPose_noz(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i)

Update pose together with VIO pose of the keyframe ignoring z axis.

Parameters
  • _T_w_i – Input translation vector3d from current pose to world.

  • _R_w_i – Input rotational matrix3d from current pose to world.

void getPoints(vector<cv::Point3f> &p_)

Get the vector of 3D landmark points of this keyframe.

Parameters

p_[out] vector of Point3f points.

void updatePoints(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i)

Update the 3D pose of all landmarks via input transform.

Parameters
  • _T_w_i – Input translational vector.

  • _R_w_i – Input rotational matrix.

void updatePoints_noz(const Eigen::Vector3d &_T_w_i, const Eigen::Matrix3d &_R_w_i)

Update the 3D pose of all landmarks via input transform, ignoring z axis.

Parameters
  • _T_w_i – Input translational vector.

  • _R_w_i – Input rotational matrix.

void reset()

Clear the loop and sequence information, only used when loading old keyframes.

void updateEnuPosition(Eigen::Vector3d &_T_w_i)

Update camera position under ENU location, only used when loading old keyframes.

Parameters

_T_w_i

void updateLoop(Eigen::Matrix<double, 8, 1> &_loop_info)

Replace loop info (relative transform) using input param.

Parameters

_loop_info

Eigen::Vector3d getLoopRelativeT()

Acquire the relative translation transform between current keyframe and its loop keyframe.

Returns

Relative translation vector3d.

double getLoopRelativeYaw()

Acquire the relative yaw angle in degree unit between current keyframe and its loop keyframe.

Returns

Yaw angle.

Eigen::Quaterniond getLoopRelativeQ()

Acquire the relative rotation quaternion between current keyframe and its loop keyframe.

Returns

Relative quaterniond.

template<class Archive>
inline void serialize(Archive &ar)

Record the variables to be serialized / de-serialized.

Template Parameters

Archive – Format of serializing (binary or XML or JSON).

Parameters

ar – The target to be serialized / de-serialized.

Public Members

double time_stamp

The keyframe creation time stamp.

int index

The keyframe unique index. For prior map case, the starting index is bigger than 1.

int local_index

Local index is only used in each time optimization. They are cleared and recalculated each time optimization is started.

Eigen::Vector3d vio_T_w_i

The current translation vector from current IMU/INS frame to initial frame.

Eigen::Matrix3d vio_R_w_i

The current rotation matrix from current IMU/INS frame to initial frame.

Eigen::Vector3d T_w_i

The current translation vector from current IMU/INS frame to world frame.

Note

Same as vio_T_w_i if no prior map is loaded. The final output is T_w_i and R_w_i.

Eigen::Matrix3d R_w_i

The current rotation matrix from current IMU/INS frame to world frame.

Note

Same as vio_T_w_i if no prior map is loaded. The final output is T_w_i and R_w_i.

Eigen::Vector3d origin_vio_T

The original VIO translation vector.

Note

If no loop detected, it is equal to vio_T_w_i.

Eigen::Matrix3d origin_vio_R

The original VIO rotation matrix.

Note

If no loop detected, it is equal to vio_R_w_i.

Eigen::Vector3d T_enu_i

The translation vector from current keyframe to ENU frame.

Note

It is only used for initial alignment. ENU frame info comes from GPS intial message.

cv::Mat image

Image of current frame for brief descriptor calculation. Released soon after that for memory efficiency.

vector<cv::Point3f> point_3d

All the 3D landmark points received from FeaturePerId::feature_per_frame output.

Note

It is calculated by feature_per

vector<cv::Point2f> point_2d_uv

2D raw points under image plane from FeaturePerId::feature_per_frame::uv output

vector<cv::Point2f> point_2d_norm

2D undistorted points under camera coordinate frame from fFeaturePerId::eature_per_frame::point output

vector<double> point_id

feature ID from FeaturePerId::feature_per_frame::feature_id output

vector<cv::KeyPoint> keypoints

Image key points in image plane generated by computeBRIEFPoint().

vector<cv::KeyPoint> keypoints_norm

Image key points in camera coordinate frame generated by computeBRIEFPoint().

vector<cv::KeyPoint> window_keypoints

Windowed key points received from point_2d_uv and generated by computeWindowBRIEFPoint().

vector<BRIEF::bitset> brief_descriptors

Key point descriptors generated by computeBRIEFPoint().

vector<BRIEF::bitset> window_brief_descriptors

Windowed key point descriptors received from point_2d_uv and generated by computeWindowBRIEFPoint().

int sequence

sequence that this keyframe belongs to (normally labeled as 1)

bool has_loop

True means this keyframe has an old keyframe loop detection.

int loop_index

If has_loop is true, loop_index means the index of that associated old keyframe.

Eigen::Matrix<double, 8, 1> loop_info

The vector containing the loop detection information.

8 elements, respectively containing 3d relative translation from this keyframe to old keyframe, 4d relative rotation quaternion, and 1d yaw angle in degree.